(!) Please ask about problems and questions regarding this tutorial on answers.ros.org. Don't forget to include in your question the link to this page, the versions of your OS & ROS, and also add appropriate tags.

Servo Controller Example

Description: Tutorial for controlling an R/C servo with rosserial and an MBED

Tutorial Level:

Next Tutorial: IR Ranger

  Show EOL distros: 

This tutorial explains how to control an R/C servo through ROS by using an MBED and rosserial. This can be used to control a release mechanism, a cheap robot arm, ROS powered biped, or anything where you need a cheap actuator. The code provided is a very basic example and shows the control of a single hobby servo.

Hardware

This example assumes that you have an MBED and a hobby r/c servo. The r/c servo can be purchased from your local hobby shop, Towerhobbies, Sparkfun, etc.

The hobby servo r/c are great little actuators because they are relatively cheap (as low as $10) but contain a gear box and motor control electronics. They are controlled by sending a squarewave pulse of 1-2 milliseconds in width every 20 milliseconds. This typically moves the servo arm from 0-180 degrees. Hobby servo's come in a huge variety of sizes, torques, and angular precision.

Code

The code for this tutorial is made extremely simple through the use of the MBED Servo library. It handles all of the low level control to generate and maintain the servo pulses. All your code needs to do is specify the pin the servo is attached to and then write the angle to the servo object. Underneath, the Servo library uses the MBED's built in timer interrupts to generate the correct pulses.

   1 /*
   2  * rosserial Servo Control Example
   3  *
   4  * This sketch demonstrates the control of hobby R/C servos
   5  * using ROS and an MBED board
   6  *
   7  */
   8 
   9 #include "mbed.h"
  10 #include "Servo.h"
  11 #include <ros.h>
  12 #include <std_msgs/UInt16.h>
  13 
  14 ros::NodeHandle  nh;
  15 
  16 #ifdef TARGET_LPC1768
  17 Servo servo(p21);
  18 #elif defined(TARGET_KL25Z) || defined(TARGET_NUCLEO_F401RE)
  19 Servo servo(D8);
  20 #else
  21 #error "You need to specify a pin for the Servo"
  22 #endif
  23 
  24 DigitalOut myled(LED1);
  25 
  26 void servo_cb( const std_msgs::UInt16& cmd_msg) {
  27     servo.position(cmd_msg.data); //set servo angle, should be from 0-180
  28     myled = !myled;  //toggle led
  29 }
  30 
  31 
  32 ros::Subscriber<std_msgs::UInt16> sub("servo", servo_cb);
  33 
  34 int main() {
  35 
  36     nh.initNode();
  37     nh.subscribe(sub);
  38 
  39     while (1) {
  40         nh.spinOnce();
  41         wait_ms(1);
  42     }
  43 }

The key servo specific areas here are the fact that we made a global Servo object, attached to the correct MBED pin, and then on every servo topic call back, we write the servos new angle to the servo object.

Testing

First, startup your roscore and the rosserial python node in their own terminal windows.

roscore

rosrun rosserial_python serial_node.py _port:=/dev/ttyACM0

rosrun rosserial_python serial_node.py /dev/ttyACM0

Now, in a new terminal window, use rostopic pub to control your servo! Simply specify the angle from 0-180 and watch it move.

rostopic pub servo std_msgs/UInt16  <angle>

Wiki: rosserial_mbed/Tutorials/Servo Controller (last edited 2015-11-20 17:22:34 by AlexisPojomovsky)